Youtube
Lie Theory 개념 정리 (SO3, SE3)
www.youtube.com
Introduction
본 포스트에서는 SLAM에서 사용되는 Lie Theory에 대해 설명한다. SLAM에서 최적화 부분을 공부하다보면 Lie Theory 기반의 최적화 방법이 자주 나오는데 해당 내용에 대한 선수지식이 없으면 최적화 과정을 이해하기 힘드므로 본 포스트에서는 SLAM의 최적화 부분을 이해하는데 필요한 핵심적인 내용을 간략하게 정리하였다. 대부분의 내용은 [6]을 참고하였다.
Group Theory
군(Group)은 집합과 두 원소의 연산인 이항 연산(binary operation)으로 이루어진 대수적 구조를 말한다. 예를 들어, 어떤 집합을
군은 일반적으로 다음과 같은 특징을 가지고 있다.
- Associativity : 군 내 임의의 세 원소
- Identity element : 군 내 임의의 원소
- Inverse : 군 내 임의의 원소
- Composition : 군 내 임의의 두 원소
Lie Group

여러 군들 중 Lie Group은 Smooth Manifold를 가지는 군을 의미한다. 이 때, Smooth Manifold란 위 그림과 같이 모든 군의 원소들이 Edge, Spike가 존재하지 않는 부드러운 상태의 Manifold를 의미하며 Lie Group은 모든 원소들이 이러한 Smooth Manifold 상에 존재하는 군을 의미한다. Smooth Manifold 상에 있는 모든 원소는 미분 가능하다는 특징이 있다.
Manifold

N차원의 Manifold
예를 들어, 임의의 quaternion

앞으로 설명할 SE(3) Lie Group의 경우는 6차원 원소가 특정 제약조건을 만족해야한다. 즉, SE(3) Lie Group의 원소는 6차원 Manifold 위에 존재해야 한다. 이는 평면 상에서 설명할 수 없으므로 3차원 구를 사용하여 설명한다.
Group Action
군의 특징 중 하나는 또 다른 집합 또는 군을 변환(=act)시킬 수 있다는 것이다. 이는 군이 특정 집합을 변환하는 연산자 역할을 할 수 있다는 것을 의미한다. 이는 Lie Theory가 3차원 공간 상에서 물체의 이동을 표현하기 적합함 도구임을 의미한다.
회전행렬
-
변환행렬
-
Topology of Lie Theory

Lie Theory의 기하학적 구조는 위 그림과 같다.
- Lie Group은 제약조건을 가지는 하나의 Manifold 상의 점들의 집합을 의미하며 non-linear한 특징을 가진다.
- Lie Algebra는 Manifold 상의 한 점인 항등원(identity element)에서 접평면(tangent space)를 의미한다. 이 때, Lie Algebra의 접평면은 오직 항등원에 접했을 때만 유효하며 linear vector space라는 특징을 가지고 있다.
Lie Group과 Lie Algebra가 중요한 이유는 두 공간 사이에 1:1 변환이 가능하기 때문이다. 따라서 복잡한 제약조건을 가진 non-linear manifold space(Lie Group)에서 연산을 직접하지 않고 비교적 간단한 linear vector space(Lie Algebra)에서 연산을 수행한 다음 이를 manifold space로 변환해주는 방식을 사용한다. 이를 가능하게 해주는 연산이 Exponential Mapping, Logarithm Mapping이다.

Exponential Mapping은 Lie Algebra → Lie Group으로 변환하는 연산을 의미하며 Logarithm Mapping은 Lie Group → Lie Algebra로 변환하는 반대의 연산을 의미한다.
Plus and Minus Operators of Lie Group
앞서 설명한 exponential mapping을 사용하면 임의의 Lie Algebra

이 때,

반대로

Tangent Space and Lie Algebra

임의의 Manifold
- 접평면
은 임의의 한 점에 대해 유일하게 결정되며 vector space이기 때문에 미적분 연산이 가능한 특징이 있다. - 접평면의 차원은 Manifold의 자유도의 개수에 의해 결정된다. 즉, SO(3)는 회전에 대한 3자유도를 가지기 때문에 so(3)는 3차원 접평면을 가지며 SE(3)는 포즈에 대한 6자유도를 가지기 때문에 se(3)는 6차원 접평면을 가진다.
- 항등원(Identity Element)에서 접평면을 특별히 Lie Algebra라고 한다.
Calculus on Lie Group

Lie Group 위에 두 원소

Jacobians on Lie Group
linear vector space에 존재하는 벡터 함수
이 때, 해당 벡터함수의 1차 편미분은 행렬이 되고 이를 특별히 자코비안(jacobian)이라고 한다.
이를 미소변화량
위와 같이 linear vector space에서는
Lie Group 상에 존재하는 벡터함수
이는 함수
자코비안

Perturbations on Lie Group
접평면이 linear vector space인 성질을 활용하여 Lie Group 원소를 확률변수의 perturbation으로 모델링 할 수 있다.

만약
이는 vector space에서 covariance의 propagataion 공식과 동일하다.
SO(3) Group

Lie Group SO(3)
SO(3) group properties
- Associativity : (
와 같이 결합 법칙이 성립한다 - Identity element :
를 만족하는 3x3 항등 행렬 이 존재한다 - Inverse :
을 만족하는 역행렬이 존재한다. 이 때 SO(3)군의 특성 상 이 된다. 즉, 이다. - Composition : SO(3)군의 합성은 아래와 같이 행렬의 곱셈 연산으로 수행한다
- Non-commutative :
교환 법칙이 성립하지 않는다 - Determinant :
을 만족한다. (Reflection, Inversion 없이 순수한 Rotation만 표현한다) - Rotation:
공간 상의 점 또는 벡터 를 다른 방향의 점 또는 벡터 로 회전시킬 수 있다. - Adjoint : 임의의 회전행렬
과 의 접평면에 존재하는 임의의 각속도 가 주어졌을 때 adjoint 행렬의 성질에 의해 다음과 같은 유용한 공식들이 도출된다.
Lie Algebra so(3)
SO(3)군의 Lie Algebra so(3)는 다음과 같은
so(3)의 생성자(Generator)들은 원점에서 각 축에 대한 회전으로부터 유도된다. 생성자는 서로 직교(orthogonal)하는 basis 행렬을 의미한다.
so(3)의 각 원소들은 생성자들의 선형결합(Linear Combination)으로 표현할 수 있다.
이 때,
Exponential Mapping and Logarithm Mapping
지수 매핑, 로그 매핑을 설명하기 앞서서 연산의 편의를 위해 일반적으로
이를 그림으로 정리하면 다음과 같다.

Lie Group SO(3)와 Lie Algebra so(3)는 지수 매핑(exponential mapping)과 로그 매핑(logarithm mapping)으로 서로 일대일 매칭되는 특징이 있다.
Exponetial Mapping의 정의에 따라
3차원 공간에서 임의의 각속도
반대칭 행렬의 특징인
가 성립한다. 위 식과 테일러 전개를 통해 식을 다시 정리하면
위 공식은 Rodrigues Formula 라고 불린다. 이는
로그 매핑은 지수 매핑의 역연산을 의미한다. 즉, 로그 매핑은 회전 행렬
-
-
만약
Derivation of Exponential Mapping
임의의 회전 행렬은 다음과 같은 성질을 만족한다.
위 식을 양측에서 시간에 대한 미분을 수행하면
이를 통해
임의의 반대칭 행렬
어떠한 반대칭 행렬에서도 그에 대응하는 벡터를 찾을 수 있다. 따라서
이 때, 방정식 왼쪽 양쪽에
시간
이 때

위 방정식은 미분방정식이므로 미분방정식의 해는 다음과 같다.
이 때,
위 식은 회전행렬이
Plus and Minus Operator of SO(3)
지금까지 설명한 exponential mapping을 사용하면 각속도

반대로

Adjoint Matrix of SO(3)

SO(3)군의 Adjoint 행렬은 임의의
각속도
so(3) 대수에 대한 Adjoint 행렬의 유도 과정은 다음과 같다.
Left and Right Jacobian of SO(3)
임의의 작은 변화량
두 방법 사이에는 다음과 같은 근사 변환 관계가 존재한다.
-
-
-
위 식에서
만약 업데이트 위치가
-
-
-
(
두 자코비안
SE(3) Group

Lie Group SE(3)
Lie 군 중 하나인 Special Euclidean 3 (SE(3))군은 3차원 공간 상에서 강체의 변환과 관련된 행렬과 이에 닫혀있는 연산들로 구성된 군을 의미한다.
SE(3) group properties
- Associativity : (
와 같이 결합 법칙이 성립한다 - Identity element :
를 만족하는 4x4 항등 행렬 이 존재한다 - Inverse :
을 만족하는 역행렬이 존재한다. - Composition : SE(3)군의 합성은 아래와 같이 행렬의 곱셈 연산으로 수행한다
- Non-commutative :
교환 법칙이 성립하지 않는다 - Transformation :
공간 상의 점 또는 벡터 를 다른 방향과 위치를 가지는 점 또는 벡터 로 변환할 수 있다.
Lie Algebra se(3)
SE(3)군의 Lie algebra se(3)는 다음과 같은
이 때,
se(3)는 다음과 같이 회전과 이동에 관련된 6개의 생성자(Generator)들이 존재한다.
se(3)의 각 원소들은 생성자들의 선형결합(Linear Combination)으로 표현할 수 있다.
Exponential Mapping and Logarithm Mapping
지수 매핑, 로그 매핑에 대해 설명하기 앞서서 SO(3)와 동일하게 연산의 편의를 위해 일반적으로
이를 그림으로 정리하면 다음과 같다.

Lie Group SE(3)와 Lie Algebra se(3)는 지수 매핑(exponential mapping)과 로그 매핑(logarithm mapping)으로 서로 일대일 매칭되는 특징이 있다. 우선, twist
se(3)의 지수 매핑은 다음과 같이 정의된다.
이 때, 회전과 관련된 부분은 SO(3)군과 동일하지만 이동과 관련된 부분은 별도의 급수 형태를 가진다.
앞서 SO(3) 파트에서 설명한 Rodrigues 공식과 반대칭 행렬의 원리를 적용하여 다시 정리하면 다음과 같다.
-
-
SE(3)군의 로그 매핑은 회전 부분은 SO(3)군의 로그 매핑을 사용하고 이동 부분은
Plus and Minus Operator of SE(3)
지금까지 설명한 exponential mapping을 사용하면 twist

반대로

Adjoint Matrix of SE(3)

SE(3)군의 Adjoint 행렬은 임의의
Twist를 다른 twist로 변환하는 행렬이므로
se(3) 대수에 대한 Adjoint 행렬의 유도 과정은 다음과 같다.
Left and Right Jacobian of SE(3)
임의의 작은 변화량
두 방법 사이에는 다음과 같은 근사 변환 관계가 존재한다.
-
-
-
-
-
위 식에서
만약 업데이트 위치가
-
-
-
-
-
(
Applications for estimation
다음으로 Lie Group을 활용한 실제 상태추정 예시를 알아본다. 아래와 같이 3차원 공간 상에 카메라와 랜드마크들이 존재한다고 가정하자.

이 때,
EKF map-based localzation

만약
카메라의 motion model과 measurement model은 다음과 같다.
-
-
이 때, 카메라의 포즈는 SE(3) 군에 속하므로
Prediction Step
-
-
Correction Step
-
위 공식은 일반적인 EKF 공식과 동일하다. 따라서 Lie Group 연산자
Pose Graph SLAM

만약
이 때, 상태변수는 다음과 같이 벡터 형태로 한 번에 묶어서 표현할 수 있다.
이 때 비선형 최적화 문제는 다음과 같이 정의할 수 있다.
이 때, residual
그리고 모든 카메라 포즈와 랜드마크에 대한 residual과 자코비안을 다음과 같이 정의할 수 있다.

위 자코비안을 활용하여 앞서 정의한 비선형 최적화 문제를 Newton step을 통해 iterative하게 풀 수 있다.
이 때 사용하는 최적화 공식 또한 Lie Group 연산자
Lie Theory-based Optimization on SLAM
3차원 공간에서 카메라 포즈를 최적화 할 때 lie group(SO(3), SE(3)) 표현법을 그대로 사용하게 되면 회전 표현법이 over-parameterized 되었기 때문에 다양한 문제점이 발생한다. over-parameterized 표현법의 단점은 다음과 같다.
- 중복되는 파라미터를 계산해야 하기 때문에 최적화 수행 시 연산량이 증가한다.
- 추가적인 자유도로 인해 수치적인 불안정성(numerical instability) 문제가 야기될 수 있다.
- 파라미터가 업데이트될 때마다 항상 제약조건을 만족하는 지 체크해줘야 한다.
반면에, lie algebra(so(3), se(3))을 사용하면 비선형 최적화(e.g., GN, LM) 방법을 통해 lie algebra의 증분량을 구하고 이를 지수 매핑 하여 lie group(SO(3), SE(3)) 공간으로 변환하면 제약조건 없는 최적화가 가능하다. 따라서 lie theory를 사용하면 기존의 constrained optimization 문제를 unconstrained opotimization 문제로 변환 하여 푸는 것과 동일한 이점이 존재한다. 또한 lie algebra는 선형 벡터공간(linear vector space)이므로 자코비안과 섭동(perturbation)을 계산하기 비교적 용이하여 기존의 최적화 기법을 적용하기 위한 모델링이 그대로 사용이 가능한 이점이 있다.

se(3) 기반 최적화를 예로 들면, SLAM에서 최적화 변수를
기존 상태의 오른쪽에 곱하느냐 왼쪽에 곱하느냐에 따라서 각각 로컬 좌표계에서 본 포즈를 업데이트할 것 인지(오른쪽) 전역 좌표계에서 본 포즈를 업데이트할 것 인지(왼쪽) 달라지게 된다.
References
1. (Paper) Lie Groups for 2D and 3D Transformations
2. (Paper) A tutorial on SE3 transformation parameterizations and on-manifold optimization
3. (Book) 입문 Visual SLAM
4. (Youtube) Modern Robotics Lecture
5. (Blog) [데이터분석] 매니폴드(manifold)란? - greatjoy
6. (Youtube) Lie theory for the roboticist (by Joan Sola)
7. (Book) State Estimation for Robotics (by Timothy Barfoot)
'Fundamental' 카테고리의 다른 글
Plücker Coordinate 개념 정리 (3) | 2022.01.05 |
---|---|
선형대수학 (Linear Algebra) 개념 정리 Part 1 (1) | 2022.01.05 |
오일러 각도 (Euler Angle) 개념 정리 (0) | 2022.01.04 |
강체 변환 (Rigid Body Transformation) 개념 정리 (0) | 2022.01.04 |
회전 행렬 (Rotation Matrix) 개념 정리 (0) | 2022.01.04 |